Skip to content


ardupilot  None  ros2  dds  micro ros  xrce  lua  sitl  scripts  plugin  gazebo  garden  SITL  debug  rangefinder  pymavlink  mavros  distance sensor  system_time  timesync  ardurover  script  cheat sheet  mavlink  wireshark  mavproxy  mission planner  cmake  gtest  ctest  101  cpp  c++  format  fmt  smart pointers  multithreading  spdlog  cyclonedds  eprosima  fastdds  aptly  apt  repository  repo  local  mirror  encryption  pgp  docker  arm  qemu  python  vscode  devcontainer  container  state  networking  network  nvidia  app  gui  tutorial  tips  volume  mount  compose  multi-stage  stage  docker compose  microsoft  dotnet  .net  c#  git  bundle  backup  submodules  github  hooks  pre-commit  marpit  presentation  marp  markdown  mermaid  mkdocs  video  ffmpeg  gstreamer  cheat-sheet  sdp  opencv  appsrc  appsink  acceleration  va-api  intel  v4l2loopback  pipe  compositor  alpha  shmsink  shmsrc  intersink  intersrc  tee  queue  udp  stream  gst  binding  gi  kml  geo  gis  spatial  gdal  ogr  raster  vector  qgc  qgroundcontrol  snippets  cheat Sheet  asyncio  event  future  thread  task  can  canbus  click  cli  cupy  numpy  gpu  dataclass  slots  dev container  fastapi  rest  uvicorn  deb  debian  package  setup  stdeb  project  jupyter  widgets  interactive  plot  matplotlib  ipywidgets  3d  subplot  open3d  point cloud  packaging  pyproject  pipx  package manager  template  black  isort  templates  cookiecutter  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  from a-z  fixture  scope  logging  pytest.ini  mock  parameterize  enum  flag  iterator  generator  yaml  yml  logging config  tuple  namedtuple  typing  annotation  generic  literal  protocol  self  typed dict  typevar  pyzmq  zmq  msgpack  slam  cartographer  slam_toolbox  build system  colcon  action  namespace  remap  control2  demo  diff-drive  ignition  ros2_control  effort  velocity  gdb  mix  multi language  qos  tag  plugins  ros  pub  sub  msg  node  time  zero-copy  shm  loan message  rmw  image  large message  discovery  zenoh  bridge  zenoh-plugin-ros2dds  algorithm  calibration  diff  pid  dev  colcon_cd  clean  custom  bloom  settings  behavior  py_trees  bt  behavior_trees  blackboard  visualization  debugging  diagnostic  DiagnosticTask  diagnostics  tutorials  math  apm  rat_runtime_monitor  bag  rosbag  rosbags  tools  smach  state machine  yasmin  web  rosbridge  vue  profile  gazebo-classic  launch  spawn  model  cook  camera  sensors  gps  imu  ray  gazebo_ros_ray_sensor  lidar  ultrsonic  range  ultrasonic  gazebo classic  wrench  gazebo_ros_state  gz  sdf  world  vscode tips  gazebogz-sim-joint-position-controller-system  simulation  ros_gz_bridge  ign  xacro  diff_drive  odom  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  tmuxp  nav  nav2  turtlebot  perception  cv_bridge  test  rclpy  goal abort  cancel goal  action client  action server  custom messages  executor  MultiThreadedExecutor  SingleThreadedExecutor  lifecycle  parameter  param  dynamic-reconfigure  get  global server  persist_parameter  service  client  setup.py  package.xml  parameters  msgs  executers  rqt  rviz  rviz2  pose  marker  tf2  local_setup  rosdep  project settings  vcstool  urdf  robot_state_publisher  urdf_to_graphiz  joint  link  robotics  path planning  trajectory  speed  filters  control  kalman_filter  kalman  filter  pcl  code  extensions  remote  ssh  json  schema  deep learning  ai  beginner  regression  reinforcement learning  q learning  gym  gymnasium  deepsort  onnx  inference  build  source  wheel  cuda  vision  siam-mask  tracking  segmentation  yolo  ultralytics  yolov8  jetson  tensorrt  rest api  js  javascript  async  cross-compiler  esp32  nano  i2c  adafruit  arduino  sensor  mb1202  uart  serial  tfmini  gpio  embedded  rpi  raspberry pi  arducam  teensy  microros  udev  rule  usb  micro python  pymakr  config  material  workshope  texture  joints  loop device  rootfs  zah  linux  rm  ubuntu  sudo  sudoers  nopasswd  visudo  shell  key  gpg  sign  commands  update-alternative  dpkg  debconf  ip  ss  netstat  snap  deploy  systemd  socat  tc  mtu  select  yocto  poky  projects  courses to follow  matrix  graphics  rotation  2d  course  drone  quad  uav  geometric control  se3  so3  joint_states  JointState  Header  vrx  buoyancy 

ROS2 update node parameter from client


Table of Content

Update parameter from other node, using set_parameters service

demo#

  • set my_int param from param basic node
terminal1: run node
ros2 run pkg_python_tutorial param_control
terminal2: list node params
ros2 param list
/basic_param:
  my_int
  use_sim_time

Know your environment#

terminal2: list node services
ros2 service list
/basic_param/describe_parameters
/basic_param/get_parameter_types
/basic_param/get_parameters
/basic_param/list_parameters
/basic_param/set_parameters
/basic_param/set_parameters_atomically
terminal2: get service interface
# get service interface
ros2 service type /basic_param/set_parameters
#
rcl_interfaces/srv/SetParameters
terminal2: show interface details
Parameter[] parameters
    string name
    ParameterValue value
        uint8 type
        bool bool_value
        int64 integer_value
        float64 double_value
        string string_value
        byte[] byte_array_value
        bool[] bool_array_value
        int64[] integer_array_value
        float64[] double_array_value
        string[] string_array_value

---
# Indicates whether setting each parameter succeeded or not and why.
SetParametersResult[] results
    bool successful
    string reason

code#

param_update_cllient.py
import rclpy
from rclpy.node import Node
from rcl_interfaces.srv import SetParameters
from rcl_interfaces.msg import Parameter, ParameterValue, ParameterType
from rcl_interfaces.srv._set_parameters import SetParameters_Response
from rcl_interfaces.msg import SetParametersResult
from rclpy.parameter_service import SetParameters

TOPIC = "/basic_param/set_parameters"

class MinimalClientAsync(Node):
    def __init__(self):
        super().__init__('update')
        self.cli = self.create_client(SetParameters, TOPIC)
        while not self.cli.wait_for_service(timeout_sec=1.0):
            self.get_logger().info('service not available, waiting again...')
        self.send_request()

    def service_call_handler(self, future):
        response: SetParameters_Response
        result: SetParametersResult
        response = future.result()
        result = response.results[0]
        self.get_logger().info(f"{result.successful}")
        self.get_logger().info(result.reason)



    def send_request(self):
        self.req = SetParameters.Request()
        param_value = ParameterValue(integer_value=150)
        param_value.type = ParameterType.PARAMETER_INTEGER
        param = Parameter(name="my_int", value=param_value)
        params = [param]
        self.req.parameters = params
        self.future = self.cli.call_async(self.req)
        self.future.add_done_callback(self.service_call_handler)

def main(args=None):
    rclpy.init(args=args)

    minimal_client = MinimalClientAsync()
    rclpy.spin(minimal_client)
    minimal_client.destroy_node()
    rclpy.shutdown()


if __name__ == "__main__":
    main()

usage#

IntRange

my_int param has limit between 10-110

terminal2
# send value 150
ros2 run pkg_python_tutorial param_update
#
[INFO] [1674974296.640533953] [update]: False
[INFO] [1674974296.640736818] [update]: Parameter my_int out of range. Min: 10, Max: 110, value: 150

# send value 100
ros2 run pkg_python_tutorial param_update
[INFO] [1674974352.207990957] [update]: True
[INFO] [1674974352.208230578] [update]

reason

set_parameters service response return SetParametersResult object for each updated parameter,
the Object has two fields
- bool successful
- string reason
When update failed reason field contain the error msg